Change MAVLink function mask back to 256 (#489)
[betaflight.git] / docs / PID tuning.md
blob932fd4277e80488d9225eff503f08af9b4795d6c
1 # PID tuning
3 Every aspect of flight dynamics is controlled by the selected "PID controller". This is an algorithm which is
4 responsible for reacting to your stick inputs and keeping the craft stable in the air by using the gyroscopes and/or
5 accelerometers (depending on your flight mode).
7 The "PIDs" are a set of tuning parameters which control the operation of the PID controller. The optimal PID settings
8 to use are different on every craft, so if you can't find someone with your exact setup who will share their settings
9 with you, some trial and error is required to find the best performing PID settings.
11 A video on how to recognise and correct different flight problems caused by PID settings is available here:
13 https://www.youtube.com/watch?v=YNzqTGEl2xQ
15 Basically, the goal of the PID controller is to bring the craft's rotation rate in all three axes to the rate that
16 you're commanding with your sticks. An error is computed which is the difference between your target rotation rate and
17 the actual one measured by the gyroscopes, and the controller tries to bring this error to zero.
19 ##PIDs
21 **The P term** controls the strength of the correction that is applied to bring the craft toward the target angle or
22 rotation rate. If the P term is too low, the craft will be difficult to control as it won't respond quickly enough to
23 keep itself stable. If it is set too high, the craft will rapidly oscillate/shake as it continually overshoots its
24 target.
26 **The I term** corrects small, long term errors. If it is set too low, the craft's attitude will slowly drift. If it is
27 set too high, the craft will oscillate (but with slower oscillations than with P being set too high).
29 **The D term** attempts to increase system stability by monitoring the rate of change in the error. If the error is rapidly converging to zero, the D term causes the strength of the correction to be backed off in order to avoid overshooting the target.
32 ##TPA and TPA Breakpoint
34 TPA stands for Throttle PID Attenuation and according to [AlexYork.net](http://blog.alexyorke.net/what-is-tpa/):
36 > "TPA basically allows an aggressively tuned multi-rotor (one that feels very locked in) to reduce its PID gains when throttle is applied beyond the TPA threshold/breakpoint in order to eliminate fast oscillations.."
38 Note that TPA is set via CLI or on the PID TUNING tab of the GUI.  tpa_breakpoint is set via CLI
40 Also note that TPA and tpa_breakpoint may not be used in certain PID Controllers.  Check the description on the individual controller.
42 TPA applies a PID value reduction in relation to full Throttle. It is used to apply dampening of PID values as full throttle is reached.
44 **TPA** = % of dampening that will occur at full throttle.
46 **tpa_breakpoint** = the point in the throttle curve at which TPA will begin to be applied.
48 An Example: With TPA = 50 (or .5 in the GUI) and tpa_breakpoint = 1500 (assumed throttle range 1000 - 2000)
50 * At 1500 on the throttle channel, the PIDs will begin to be dampened.
51 * At 3/4 throttle (1750), PIDs are reduced by approximately 25% (half way between 1500 and 2000 the dampening will be 50% of the total TPA value of 50% in this example)
52 * At full throttle (2000) the full amount of dampening set in TPA is applied. (50% reduction in this example)
53 * TPA can lead into increase of rotation rate when more throttle applied. You can get faster flips and rolls when more throttle applied due to coupling of PID's and rates. Only PID controllers MWREWRITE and LUX are using linear TPA implementation, where no rotation rates are affected when TPA is being used.
55 ![tpa example chart](https://cloud.githubusercontent.com/assets/1668170/6053290/655255dc-ac92-11e4-9491-1a58d868c131.png "TPA Example Chart")
58 **How and Why to use this?**
60 If you are getting oscillations starting at say 3/4 throttle, set tpa breakpoint = 1750 or lower (remember, this is assuming your throttle range is 1000-2000), and then slowly increase TPA until your oscillations are gone. Usually, you will want tpa breakpoint to start a little sooner then when your oscillations start so you'll want to experiment with the values to reduce/remove the oscillations.
62 ## PID controllers
64 INAV has 3 built-in PID controllers which each have different flight behavior. Each controller requires
65 different PID settings for best performance, so if you tune your craft using one PID controller, those settings will
66 likely not work well on any of the other controllers.
68 You can change between PID controllers by running `set pid_controller=x` on the CLI tab of the INAV
69 Configurator, where `x` is the controller you want to use. Please read these notes first before trying one
70 out.
72 Note that older INAV versions had 6 pid controllers, experimental and old ones were removed in 1.11.0 / API 1.14.0.
74 ### PID controller "MW23"
76 This PID Controller is a direct port of the PID controller from MultiWii 2.3 and later.
78 The algorithm is handling roll and pitch differently to yaw. Users with problems on yaw authority should try this one.
80 In Horizon and Angle modes, this controller uses both the LEVEL "P" and "I" settings in order to tune the
81 auto-leveling corrections in a similar way to the way that P and I settings are applied to roll and yaw axes in the acro
82 flight modes. The LEVEL "D" term is used as a limiter to constrain the maximum correction applied by the LEVEL "P" term.
84 ### PID controller "MWREWRITE"
86 This is a newer PID controller that is derived from the one in MultiWii 2.3 and later. It works better from
87 all accounts, and fixes some inherent problems in the way the old one worked. From reports, tuning is apparently easier,
88 and it tolerates a wider range of PID values well.
90 In Angle mode, this controller uses the LEVEL "P" PID setting to decide how strong the auto-level correction should
91 be. Note that the default value for P_Level is 90.  This is more than likely too high of a value for most, and will cause the model to be very unstable in Angle Mode, and could result in loss of control.  It is recommended to change this value to 20 before using PID Controller 1 in Angle Mode.
93 In Horizon mode, this controller uses the LEVEL "I" PID setting to decide how much auto-level correction should be applied. Level "I" term: Strength of horizon auto-level. value of 0.030 in the configurator equals to 3.0 for Level P. Level "D" term: Strength of horizon transition. 0 is more stick travel on level and 255 is more rate mode what means very narrow angle of leveling.
95 ### PID controller "LUX"
97 This is a new floating point based PID controller. MW23 and MWREWRITE use integer arithmetic, which was faster in the days of the
98 slower 8-bit MultiWii controllers, but is less precise.
100 This controller has code that attempts to compensate for variations in the looptime, which should mean that the PIDs
101 don't have to be retuned when the looptime setting changes.
103 There were initially some problems with horizon mode, and sluggishness in acro mode, that were recently fixed by
104 nebbian in v1.6.0.
106 It is the first PID Controller designed for 32-bit processors and not derived from MultiWii.
108 The strength of the auto-leveling correction applied during Angle mode is set by the parameter "level_angle" which
109 is labeled "LEVEL Proportional" in the GUI. This can be used to tune the auto-leveling strength in Angle mode compared to
110 Horizon mode. The default is 5.0.
112 The strength of the auto-leveling correction applied during Horizon mode is set by the parameter "level_horizon" which
113 is labeled "LEVEL Integral" in the GUI. The default is 3.0, which makes the Horizon mode apply weaker self-leveling than
114 the Angle mode. Note: There is currently a bug in the Configurator which shows this parameter divided by 100 (so it
115 shows as 0.03 rather than 3.0).
117 The transition between self-leveling and acro behavior in Horizon mode is controlled by the "sensitivity_horizon"
118 parameter which is labeled "LEVEL Derivative" in the INAV Configurator GUI. This sets the percentage of your
119 stick travel that should have self-leveling applied to it, so smaller values cause more of the stick area to fly using
120 only the gyros. The default is 75%
122 For example, at a setting of "100" for "sensitivity_horizon", 100% self-leveling strength will be applied at center
123 stick, 50% self-leveling will be applied at 50% stick, and no self-leveling will be applied at 100% stick. If
124 sensitivity is decreased to 75, 100% self-leveling will be applied at center stick, 50% will be applied at 63%
125 stick, and no self-leveling will be applied at 75% stick and onwards.
127 ## RC rate, Pitch and Roll Rates (P/R rate before they were separated), and Yaw rate
129 ### RC Rate
131 An overall multiplier on the RC stick inputs for pitch, rol;, and yaw.
133 On PID Controller MW23 can be used to set the "feel" around center stick for small control movements. (RC Expo also affects this).For PID Controllers MWREWRITE and LUX, this basically sets the baseline stick sensitivity
135 ### Pitch and Roll rates
137 In PID Controller MW23 the affect of the PID error terms for P and D are gradually lessened as the control sticks are moved away from center, ie 0.3 rate gives a 30% reduction of those terms at full throw, effectively making the stabilizing effect of the PID controller less at stick extremes. This results in faster rotation rates. So for these controllers, you can set center stick sensitivity to control movement with RC rate above, and yet have much faster rotation rates at stick extremes.
139 For PID Controllers MWREWRITE and LUX, this is an multiplier on overall stick sensitivity, like RC rate, but for roll and pitch independently. Stablility (to outside factors like turbulence) is not reduced at stick extremes. A zero value is no increase in stick sensitivity over that set by RC rate above. Higher values increases stick sensitivity across the entire stick movement range.
141 ### Yaw Rate
143 In PID Controllers MWREWRITE and LUX, it acts as a stick sensitivity multiplier, as explained above.